Using a ROS Node

You can update the controller parameters from your node. Here is a simple example:

   1 import roslib; roslib.load_manifest('sr_hand')
   2 import rospy
   3 
   4 from sr_robot_msgs.msg import joint, sendupdate, contrlr
   5 
   6 def talker():
   7     pub2 = rospy.Publisher('contrlr', contrlr)
   8     data_to_send = ["p:0","i:0"]
   9     pub2.publish( contrlr( contrlr_name="smart_motor_ff2" , 
  10                            list_of_parameters = data_to_send, 
  11                            length_of_list = len(data_to_send) ) )
  12 
  13 if __name__ == '__main__':
  14     try:
  15         talker()
  16     except rospy.ROSInterruptException: pass

In the data_to_send vector, you have a list of possible parameters you can modify. The description of those parameters is made in the standard doc you received with the hardware, describing them is out of the scope for this tutorial.

  • int16 p
  • int16 i
  • int16 d
  • int16 imax
  • int16 target
  • int16 sensor
  • int16 valve
  • int16 deadband
  • int16 offset
  • int16 shift
  • int16 max
  • int16 motor_maxforce
  • int16 motor_safeforce
  • int16 force_p
  • int16 force_i
  • int16 force_d
  • int16 force_imax
  • int16 force_out_shift
  • int16 force_deadband
  • int16 force_offset
  • int16 sensor_imax
  • int16 sensor_deadband
  • int16 sensor_offset
  • int16 max_temperature
  • int16 max_current

Using the Command Line

You can publish the contrlr message using rostopic:

$ rostopic pub /srh/contrlr sr_robot_msgs/contrlr "{contrlr_name: smart_motor_ff2, list_of_parameters: [\"p:0\",\"i:0\"], length_of_list: 1}"

Wiki: sr_hand/Tutorialcontent/Setting new Controller Parameters Electric (last edited 2013-05-03 07:01:07 by AndrewPether)